Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags. |
Train objects from bagfiles
Description: Learn how to train object models form bagfiles given by the 'solution in perception challenge' datasetKeywords: object training, Care-O-bot
Tutorial Level: INTERMEDIATE
Train from bagfiles
Record Image Process
Run cob_object_detection
roslaunch cob_object_detection object_detection.launch
cob_object_detection will assume the presence of the following topics within the bagfiles
color image <sensor_msgs::Image>
point cloud <sensor_msgs::PointCloud2>
object pose <cob_object_detection_msgs::PoseRT>
color image mask <sensor_msgs::Image>
camera info <sensor_msgs::CameraInfo>
Before you play the bagfile you have to assign an object name to the dataset, either by using dynamic reconfigure
rosrun dynamic_reconfigure reconfigure_gui
or by using a ROS servicecall
rosservice call /object_detection/train_object_rename_bagfile ["obj_01"]
Now, you are ready to play the bagfiles, with "-r" option to lower the speed in order to prevent topics from being dropped.
rosbag play <file> -r 0.3
cob_object_detection synchronises the images and converts the training data to the cob_object_detection specific file format.
Build models
After recording the data you can build an object model by calling
rosservice call /object_detection/train_object_bagfile ["<object name>"]
Detect from bagfiles
In order to test the detection of the trained models on the bagfiles, launch cob_object_detection (if not already running) and make that all objects are loaded.
roslaunch cob_object_detection object_detection.launch
Then play the bagfile.
rosbag play <file>
cob_object_detection will synchronise with the topics:
color image <sensor_msgs::Image>
point cloud <sensor_msgs::PointCloud2>
pose <geometry_msgs::PoseStamped>
Camera Info <sensor_msgs::CameraInfo>
You can compare the detection results with the object mapping from the bagefile. Each Object is positioned in a predefined slot.
Test Data
Test data is available at solution in perception challenge website, or directly here